Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

AP_Relay: Refactor to support RELAYx_FUNCTION #25108

Merged
merged 16 commits into from
Dec 18, 2023

Conversation

WickedShell
Copy link
Contributor

@WickedShell WickedShell commented Sep 26, 2023

This refactors the AP_Relay library as proposed on the dev call yesterday.

Things that stand out from the refactoring:

  • You can now have per pin defaults. This is something I've been desperate for, because a number of our devices need opposite polarity. I've actually handled this in the past with inverters, but it's still frustrating.
  • Each relay is hidden as an enable parameter, so you don't see/notice the cost of the extra default/function parameters unless you are using a given relay
  • There was a small edge case before where changing a pair of relays one after the other (such as what we have to do in ICE), would result in logging just the first change, this now will catch both of these, but still rate limits logging.
  • In order to walk through the parameters, you need to have an update call, but this is part of what made the logging handling above better.
  • If a relay has a key feature assigned to it (say in this case ignition), a GCS user can't accidentally send the wrong relay command and turn off their ignition. This is actually a very significant win for my use cases. I have some relay outputs that scripts currently control, and the user has been known to try and toggle them with the relay interface in MP, which has resulted in very erroneous (and semi dangerous output). If we add some scripting functions to the list this entire failure mode disappears.

Downsides:

  • If you are using all 6 relays then you will be viewing more parameters then before. As we start to refactor away various libraries to use this interface we should see that reduced.
  • Initial setup is a bit more complicated because changing the function is an enable parameter, necessitating a param download.

Things missing as currently presented:

  • Parameter conversion
  • Need to correct that the params currently show up as RELAY_X_FUNCTION and the like. That's straightforward.

I haven't done the work to do parameter conversion yet, I wanted to present a prototype that is working with a CubeOrangePlus on the bench, with a oscilloscope hooked up to the outputs. Pin states were toggled using both the relay and engine commands in MAVProxy.

@magicrub magicrub changed the title AP_Relay: Refactor to support RELAYX_FUNCTION AP_Relay: Refactor to support RELAYx_FUNCTION Sep 26, 2023
@Hwurzburg Hwurzburg added the WikiNeeded needs wiki update label Sep 27, 2023
libraries/AP_Relay/AP_Relay_Params.cpp Outdated Show resolved Hide resolved
@WickedShell WickedShell marked this pull request as ready for review October 4, 2023 00:18
libraries/AP_Relay/AP_Relay_Params.cpp Outdated Show resolved Hide resolved
// @User: Standard
AP_GROUPINFO("PIN", 2, AP_Relay_Params, pin, -1),

// @Param: DEFAULT
Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

what is the state during boot period for a pin that will become a relay output?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It's defined by the hwdef (both bootloader and normal firmware) + any hardware level pullups. This is the same as it always has been, and there is no provision to let you control the pins from the bootloader.

tridge
tridge previously requested changes Oct 23, 2023
Copy link
Contributor

@tridge tridge left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we should try to remove the update() call, and do the logging at the time the set or toggle, to avoid excessive logging we will need a hal.gpio read first so we only log when the value actually changes
also removing _pin_states will avoid race conditions

libraries/AP_Relay/AP_Relay_Params.h Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.h Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
@WickedShell
Copy link
Contributor Author

I think we should try to remove the update() call, and do the logging at the time the set or toggle, to avoid excessive logging we will need a hal.gpio read first so we only log when the value actually changes
also removing _pin_states will avoid race conditions

Done. Generally it's more readable (although with comments it didn't end up shorter). The only thing I'm aware of is that when you start logging you might not get any indication of where a relay was before you started. And sending out the MAVLink message requires scanning all the pins.

@tridge
Copy link
Contributor

tridge commented Nov 13, 2023

@WickedShell we can't really do anything on the dev call with it failing the relay CI tests. Did you want someone else to work on it?

@rmackay9
Copy link
Contributor

looking forward to this restructure.

Copy link
Contributor

@rmackay9 rmackay9 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

Copy link
Contributor

@peterbarker peterbarker left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Looks fine, really.

Has the Rover change been tested in SITL?

Tools/autotest/rover.py Outdated Show resolved Hide resolved
} else {
ap_relay->on(0);
}
ap_relay->set(AP_Relay_Params::FUNCTION::CAMERA, !_params.relay_on);
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This pattern precludes us having two relay cameras, it seems. You might be in the second camera backend here.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Your right, but this is the current behavior. We certainly could add a second camera relay function in the future.

libraries/AP_Parachute/AP_Parachute.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay.cpp Outdated Show resolved Hide resolved
libraries/AP_Relay/AP_Relay_Params.h Outdated Show resolved Hide resolved
Tools/autotest/arduplane.py Outdated Show resolved Hide resolved
@IamPete1
Copy link
Member

Has the Rover change been tested in SITL?

Yes, tested param conversion and arming check in SITL. I have not tested the actual relay outputs, but CI covers lots of the other functions.

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

7 participants